Skip to content


ai  101  pytorch  classification  nvidia  cuda  install  tensorrt  yolo  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  cmake  gtest  ctest  cpp  c++  format  fmt  multithreading  spdlog  camera  coordinate system  orb  matching  opencv  build  transformation  computer vision  homography  optical flow  of  trackers  cv  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  tips  ign-transport  sensors  lidar  aptly  apt  encryption  pgp  docker  git  bundle  github  hooks  pre-commit  lxd  container  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  snippets  cheat Sheet  python  asyncio  future  click  cli  numpy  project  template  black  isort  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  mock  iterator  generator  logging  tuple  namedtuple  typing  annotation  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  gdb  qos  tag  plugins  msg  node  zero-copy  shm  tutorial  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  rpi  arm  qemu  settings  behavior  plot  visualization  debugging  diagnostic  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  effort  odom  ign  gz  xacro  ros_ign  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  deb  package  setup  local_setup  rosdep  package manager  project settings  vcstool  cross-compiler  nano  texture  tmuxp  rootfs  embedded  zah  linux  rm  ubuntu  udev  ip  ss  network  netstat  snap  deploy  ssh  systemd  mkdocs  extensions  socat  networking  serial  udp  tc  mtu  select  px4  robotics  kalman_filter  kalman  filter  control  todo  vscode-ext  json  yaml  schema  yocto  poky  world  gazebo_ros2_control  position_controller  effort_controller  velocity_controller  urdf  gazebo_ros_force  gazebo_ros_joint_state_publisher  robot_state_publisher  joint_state_publisher  projects  vrx  buoyancy 

ROS2 update node parameter from client


Table of Content

Update parameter from other node, using set_parameters service

demo#

  • set my_int param from param basic node
terminal1: run node
ros2 run pkg_python_tutorial param_control
terminal2: list node params
ros2 param list
/basic_param:
  my_int
  use_sim_time

Know your environment#

terminal2: list node services
ros2 service list
/basic_param/describe_parameters
/basic_param/get_parameter_types
/basic_param/get_parameters
/basic_param/list_parameters
/basic_param/set_parameters
/basic_param/set_parameters_atomically
terminal2: get service interface
# get service interface
ros2 service type /basic_param/set_parameters
#
rcl_interfaces/srv/SetParameters
terminal2: show interface details
Parameter[] parameters
    string name
    ParameterValue value
        uint8 type
        bool bool_value
        int64 integer_value
        float64 double_value
        string string_value
        byte[] byte_array_value
        bool[] bool_array_value
        int64[] integer_array_value
        float64[] double_array_value
        string[] string_array_value

---
# Indicates whether setting each parameter succeeded or not and why.
SetParametersResult[] results
    bool successful
    string reason

code#

param_update_cllient.py
import rclpy
from rclpy.node import Node
from rcl_interfaces.srv import SetParameters
from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType
from rcl_interfaces.srv._set_parameters import SetParameters_Response
from rcl_interfaces.msg import SetParametersResult
from rclpy.parameter_service import SetParameters

TOPIC = "/basic_param/set_parameters"

class MinimalClientAsync(Node):
    def __init__(self):
        super().__init__('update')
        self.cli = self.create_client(SetParameters, TOPIC)
        while not self.cli.wait_for_service(timeout_sec=1.0):
            self.get_logger().info('service not available, waiting again...')
        self.send_request()

    def service_call_handler(self, future):
        response: SetParameters_Response
        result: SetParametersResult
        response = future.result()
        result = response.results[0]
        self.get_logger().info(f"{result.successful}")
        self.get_logger().info(result.reason)



    def send_request(self):
        self.req = SetParameters.Request()
        param_value = ParameterValue(integer_value=150)
        param_value.type = ParameterType.PARAMETER_INTEGER
        param = Parameter(name="my_int", value=param_value)
        params = [param]
        self.req.parameters = params
        self.future = self.cli.call_async(self.req)
        self.future.add_done_callback(self.service_call_handler)

def main(args=None):
    rclpy.init(args=args)

    minimal_client = MinimalClientAsync()
    rclpy.spin(minimal_client)
    minimal_client.destroy_node()
    rclpy.shutdown()


if __name__ == "__main__":
    main()

usage#

IntRange

my_int param has limit between 10-110

terminal2
# send value 150
ros2 run pkg_python_tutorial param_update
#
[INFO] [1674974296.640533953] [update]: False
[INFO] [1674974296.640736818] [update]: Parameter my_int out of range. Min: 10, Max: 110, value: 150

# send value 100
ros2 run pkg_python_tutorial param_update
[INFO] [1674974352.207990957] [update]: True
[INFO] [1674974352.208230578] [update]

reason

set_parameters service response return SetParametersResult object for each updated parameter,
the Object has two fields
- bool successful
- string reason
When update failed reason field contain the error msg